Skip to content

Conversation

@sloretz
Copy link
Contributor

@sloretz sloretz commented Jul 25, 2022

This enables the TFListener to get the authority, that is the name of the node containing the publisher who published the transform.

This doesn't enable tf2_monitor to get the authority. I didn't see a good API to get the data there, so I left it unresolved.

@sloretz sloretz added the enhancement New feature or request label Jul 25, 2022
@sloretz sloretz self-assigned this Jul 25, 2022
@sloretz
Copy link
Contributor Author

sloretz commented Jul 25, 2022

CI (build: --packages-above-and-dependencies tf2_ros test: --packages-above tf2_ros)

  • Linux Build Status
  • Linux-aarch64 Build Status
  • Windows Build Status


TEST(transform_listener, authority_present)
{
const std::string pub_namespace = "/tflistnertest/ns";
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
const std::string pub_namespace = "/tflistnertest/ns";
const std::string pub_namespace = "/tflistenertest/ns";

auto listener = tf2_ros::TransformListener(buffer, listener_node);

// Wait for pub/sub to match
while(pub->get_subscription_count() == 0) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
while(pub->get_subscription_count() == 0) {
while (pub->get_subscription_count() == 0) {

Also, can we put a timeout on this? In case this fails for some reason, I'd prefer this didn't hang forever.

pub->publish(msg);

// Wait for sub to get message
while(!buffer.canTransform("parent", "child", tf2::TimePointZero)) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Suggested change
while(!buffer.canTransform("parent", "child", tf2::TimePointZero)) {
while (!buffer.canTransform("parent", "child", tf2::TimePointZero)) {

Same comment here about adding a timeout.

Comment on lines +82 to +84
const std::string as_yaml = buffer.allFramesAsYAML();
EXPECT_TRUE(as_yaml.find(pub_node_name) != std::string::npos) << as_yaml;
EXPECT_TRUE(as_yaml.find(pub_namespace) != std::string::npos) << as_yaml;
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I know that this is the easiest way to do this, but it seems imprecise. That is, we aren't really checking that the authority was set properly; we're just checking whether the node name exists anywhere in that YAML, which could happen for other reasons. Is there a way we could make these checks more precise?

Comment on lines +77 to +80
for (const rclcpp::TopicEndpointInfo & pub : endpoints) {
// Compare gid to see if this is the right publisher
bool match = true;
for (decltype(RMW_GID_STORAGE_SIZE) i = 0; i < RMW_GID_STORAGE_SIZE; ++i) {
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'm somewhat concerned about the performance impact of this check, particularly on networks with lots of /tf publishers. While I know that the inner loop has a fixed number of iterations, it is still the case that we are going to be doing this linear search on every single reception of a tf2 frame, which seems expensive. Should we consider a map or an unordered_map here?

Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

@clalancette you mean, keeping an updated map GID -> EndpointInfo, in order to simplify this part of code by retrieving the node by key GID?

std::unordered_map would be a good choice? What are the numerical properties of Node GIDs? Are there known specific/custom hashing strategies used somewhere else to take into account?

I'm trying to figure out what this one needs to get merged. Other comments seem easy fixes.

_make_authority_str(
const std::vector<rclcpp::TopicEndpointInfo> & endpoints,
const rmw_gid_t & pub_gid,
std::string & authority)
Copy link
Contributor

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is a nit, but instead of an output authority variable, maybe we can have this function return std::string, with an empty string meaning "not found"? I'm not sure if that API is better, so feel free to disregard this comment if you don't like it.

@clalancette
Copy link
Contributor

@sloretz What is the status of this PR? Do you think you might pick it back up, or should we close it for now?

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

enhancement New feature or request

Projects

None yet

Development

Successfully merging this pull request may close these issues.

4 participants